From 98ba554fdcf1b59d3f948fb673391ee6b0162847 Mon Sep 17 00:00:00 2001 From: Shingo Matsuura Date: Sun, 6 Nov 2016 09:42:19 +0900 Subject: [PATCH] AP_RangeFinder: change comment about fall through LEDDARONE_MODBUS_INIT case --- libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index 37c9d7fd78..483ac126ee 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -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