From 1ffd69776915daa3fc6a2ff642118570a8c7e7c0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Jan 2020 20:12:06 +1100 Subject: [PATCH] Copter: add missing fallthrough statements --- ArduCopter/mode_althold.cpp | 2 +- ArduCopter/mode_flowhold.cpp | 2 +- ArduCopter/mode_loiter.cpp | 2 +- ArduCopter/mode_poshold.cpp | 2 +- ArduCopter/mode_sport.cpp | 2 +- ArduCopter/mode_stabilize_heli.cpp | 1 + 6 files changed, 6 insertions(+), 5 deletions(-) diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 548a918c41..ecd0b5d1b9 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -55,7 +55,7 @@ void ModeAltHold::run() case AltHold_Landed_Ground_Idle: attitude_control->set_yaw_target_to_current_heading(); - // FALLTHROUGH + FALLTHROUGH; case AltHold_Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms(); diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index ab92a8242b..1bd4e244e1 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -283,7 +283,7 @@ void ModeFlowHold::run() case AltHold_Landed_Ground_Idle: attitude_control->set_yaw_target_to_current_heading(); - // FALLTHROUGH + FALLTHROUGH; case AltHold_Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms(); diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 8597624c14..b62233513e 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -151,7 +151,7 @@ void ModeLoiter::run() case AltHold_Landed_Ground_Idle: attitude_control->set_yaw_target_to_current_heading(); - // FALLTHROUGH + FALLTHROUGH; case AltHold_Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms(); diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index cc4e435e91..676d3faea3 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -150,7 +150,7 @@ void ModePosHold::run() loiter_nav->init_target(); loiter_nav->update(); attitude_control->set_yaw_target_to_current_heading(); - // FALLTHROUGH + FALLTHROUGH; case AltHold_Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms(); diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 0b0fa1f51d..f411424b67 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -103,7 +103,7 @@ void ModeSport::run() case AltHold_Landed_Ground_Idle: attitude_control->set_yaw_target_to_current_heading(); - // FALLTHROUGH + FALLTHROUGH; case AltHold_Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms(); diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index 633d0396c0..93029ea346 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -65,6 +65,7 @@ void ModeStabilize_Heli::run() if (!motors->limit.throttle_lower) { set_land_complete(false); } + break; case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::SPOOLING_DOWN: // do nothing