Browse Source

AP_Radio: fix fallthrough with ArduPilot macro

master
Pierre Kancir 7 years ago committed by Francisco Ferreira
parent
commit
43c6f87290
  1. 2
      libraries/AP_Radio/AP_Radio_cc2500.cpp
  2. 4
      libraries/AP_Radio/AP_Radio_cypress.cpp

2
libraries/AP_Radio/AP_Radio_cc2500.cpp

@ -573,7 +573,7 @@ void AP_Radio_cc2500::irq_handler(void) @@ -573,7 +573,7 @@ void AP_Radio_cc2500::irq_handler(void)
case STATE_SEARCH:
protocolState = STATE_DATA;
// fallthrough
FALLTHROUGH;
case STATE_DATA: {
bool ok = false;

4
libraries/AP_Radio/AP_Radio_cypress.cpp

@ -1138,7 +1138,7 @@ void AP_Radio_cypress::irq_handler(void) @@ -1138,7 +1138,7 @@ void AP_Radio_cypress::irq_handler(void)
switch (state) {
case STATE_AUTOBIND:
// fallthrough
FALLTHROUGH;
case STATE_RECV:
case STATE_BIND:
irq_handler_recv(rx_status);
@ -1191,7 +1191,7 @@ void AP_Radio_cypress::irq_timeout(void) @@ -1191,7 +1191,7 @@ void AP_Radio_cypress::irq_timeout(void)
case STATE_AUTOBIND:
case STATE_SEND_TELEM_WAIT:
state = STATE_RECV;
// fall through
FALLTHROUGH;
default:
write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END);
write_register(CYRF_RX_ABORT, 0);

Loading…
Cancel
Save