Copter: add missing fallthrough statements

This commit is contained in:
Peter Barker 2020-01-09 20:12:06 +11:00 committed by Peter Barker
parent f6bb94ff33
commit 1ffd697769
6 changed files with 6 additions and 5 deletions

View File

@ -55,7 +55,7 @@ void ModeAltHold::run()
case AltHold_Landed_Ground_Idle: case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH FALLTHROUGH;
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();

View File

@ -283,7 +283,7 @@ void ModeFlowHold::run()
case AltHold_Landed_Ground_Idle: case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH FALLTHROUGH;
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();

View File

@ -151,7 +151,7 @@ void ModeLoiter::run()
case AltHold_Landed_Ground_Idle: case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH FALLTHROUGH;
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();

View File

@ -150,7 +150,7 @@ void ModePosHold::run()
loiter_nav->init_target(); loiter_nav->init_target();
loiter_nav->update(); loiter_nav->update();
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH FALLTHROUGH;
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();

View File

@ -103,7 +103,7 @@ void ModeSport::run()
case AltHold_Landed_Ground_Idle: case AltHold_Landed_Ground_Idle:
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
// FALLTHROUGH FALLTHROUGH;
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();

View File

@ -65,6 +65,7 @@ void ModeStabilize_Heli::run()
if (!motors->limit.throttle_lower) { if (!motors->limit.throttle_lower) {
set_land_complete(false); set_land_complete(false);
} }
break;
case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN: case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing // do nothing