Browse Source

Copter: add missing fallthrough statements

c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
1ffd697769
  1. 2
      ArduCopter/mode_althold.cpp
  2. 2
      ArduCopter/mode_flowhold.cpp
  3. 2
      ArduCopter/mode_loiter.cpp
  4. 2
      ArduCopter/mode_poshold.cpp
  5. 2
      ArduCopter/mode_sport.cpp
  6. 1
      ArduCopter/mode_stabilize_heli.cpp

2
ArduCopter/mode_althold.cpp

@ -55,7 +55,7 @@ void ModeAltHold::run() @@ -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();

2
ArduCopter/mode_flowhold.cpp

@ -283,7 +283,7 @@ void ModeFlowHold::run() @@ -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();

2
ArduCopter/mode_loiter.cpp

@ -151,7 +151,7 @@ void ModeLoiter::run() @@ -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();

2
ArduCopter/mode_poshold.cpp

@ -150,7 +150,7 @@ void ModePosHold::run() @@ -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();

2
ArduCopter/mode_sport.cpp

@ -103,7 +103,7 @@ void ModeSport::run() @@ -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();

1
ArduCopter/mode_stabilize_heli.cpp

@ -65,6 +65,7 @@ void ModeStabilize_Heli::run() @@ -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

Loading…
Cancel
Save