mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 09:53:58 -04:00
AP_RangeFinder: use FALLTHROUGH define
When falling through on a case switch, allow to add an empty statement with the correct attribute to tell the compiler this behavior is intended.
This commit is contained in:
parent
b37ca322f1
commit
7b0d6166e1
@ -71,14 +71,17 @@ bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
|
|||||||
read_len = 0;
|
read_len = 0;
|
||||||
modbus_status = LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST;
|
modbus_status = LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST;
|
||||||
}
|
}
|
||||||
// no break to fall through to next state LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST immediately
|
|
||||||
|
// fall through to next state LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST
|
||||||
|
// immediately
|
||||||
|
FALLTHROUGH;
|
||||||
|
|
||||||
case LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST:
|
case LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST:
|
||||||
// send a request message for Modbus function 4
|
// send a request message for Modbus function 4
|
||||||
uart->write(send_request_buffer, sizeof(send_request_buffer));
|
uart->write(send_request_buffer, sizeof(send_request_buffer));
|
||||||
modbus_status = LEDDARONE_MODBUS_STATE_SENT_REQUEST;
|
modbus_status = LEDDARONE_MODBUS_STATE_SENT_REQUEST;
|
||||||
last_sending_request_ms = AP_HAL::millis();
|
last_sending_request_ms = AP_HAL::millis();
|
||||||
// no break
|
FALLTHROUGH;
|
||||||
|
|
||||||
case LEDDARONE_MODBUS_STATE_SENT_REQUEST:
|
case LEDDARONE_MODBUS_STATE_SENT_REQUEST:
|
||||||
if (uart->available()) {
|
if (uart->available()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user