mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: add missing fallthrough statements
This commit is contained in:
parent
f6bb94ff33
commit
1ffd697769
@ -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();
|
||||||
|
@ -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();
|
||||||
|
@ -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();
|
||||||
|
@ -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();
|
||||||
|
@ -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();
|
||||||
|
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user