diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index cd191397404ebd..2af836a45542fc 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -56,16 +56,14 @@ void ModeAcro_Heli::run() attitude_control->reset_rate_controller_I_terms_smoothly(); } break; + case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + case AP_Motors::SpoolState::SPOOLING_DOWN: if (copter.ap.land_complete && !motors->using_leaky_integrator()) { attitude_control->reset_target_and_rate(false); attitude_control->reset_rate_controller_I_terms_smoothly(); } break; - case AP_Motors::SpoolState::SPOOLING_UP: - case AP_Motors::SpoolState::SPOOLING_DOWN: - // do nothing - break; } if (!motors->has_flybar()){ diff --git a/ArduCopter/mode_drift.cpp b/ArduCopter/mode_drift.cpp index 2897015f03b2df..3cf53551f86ca3 100644 --- a/ArduCopter/mode_drift.cpp +++ b/ArduCopter/mode_drift.cpp @@ -106,7 +106,9 @@ void ModeDrift::run() } break; + case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + case AP_Motors::SpoolState::SPOOLING_DOWN: // clear landing flag above zero throttle if (!copter.is_tradheli()) { if (!motors->limit.throttle_lower) { @@ -119,11 +121,6 @@ void ModeDrift::run() } } break; - - case AP_Motors::SpoolState::SPOOLING_UP: - case AP_Motors::SpoolState::SPOOLING_DOWN: - // do nothing - break; } // call attitude controller diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index 00cf7eb47df158..20dccc5b964b30 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -63,16 +63,14 @@ void ModeStabilize_Heli::run() attitude_control->reset_rate_controller_I_terms_smoothly(); } break; + case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + case AP_Motors::SpoolState::SPOOLING_DOWN: if (copter.ap.land_complete && !motors->using_leaky_integrator()) { attitude_control->reset_target_and_rate(false); attitude_control->reset_rate_controller_I_terms_smoothly(); } break; - case AP_Motors::SpoolState::SPOOLING_UP: - case AP_Motors::SpoolState::SPOOLING_DOWN: - // do nothing - break; } // call attitude controller