diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 3af360a1df..732e8f1a8f 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -27,7 +27,7 @@ void ModeAcro::run() switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: // Motors Stopped - attitude_control->reset_target_and_rate(); + attitude_control->reset_target_and_rate(true); attitude_control->reset_rate_controller_I_terms(); break; diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index 89f256c2f6..6c9a2b967c 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -45,14 +45,14 @@ void ModeAcro_Heli::run() switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: // Motors Stopped - attitude_control->reset_target_and_rate(); + attitude_control->reset_target_and_rate(false); attitude_control->reset_rate_controller_I_terms(); break; case AP_Motors::SpoolState::GROUND_IDLE: // If aircraft is landed, set target heading to current and reset the integrator // Otherwise motors could be at ground idle for practice autorotation if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) { - attitude_control->reset_target_and_rate(); + attitude_control->reset_target_and_rate(false); attitude_control->reset_rate_controller_I_terms_smoothly(); } break; diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index b272cdd823..a1e303f485 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -50,7 +50,7 @@ void ModeAltHold::run() case AltHold_MotorStopped: attitude_control->reset_rate_controller_I_terms(); - attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; diff --git a/ArduCopter/mode_drift.cpp b/ArduCopter/mode_drift.cpp index 752727cf9a..bfd85ed4be 100644 --- a/ArduCopter/mode_drift.cpp +++ b/ArduCopter/mode_drift.cpp @@ -91,7 +91,7 @@ void ModeDrift::run() switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: // Motors Stopped - attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_yaw_target_and_rate(false); attitude_control->reset_rate_controller_I_terms(); break; diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index d43dfb386a..b6e031bf66 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -102,7 +102,7 @@ void ModePosHold::run() case AltHold_MotorStopped: attitude_control->reset_rate_controller_I_terms(); - attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 9051c97eb8..1763c3df33 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -76,7 +76,7 @@ void ModeSport::run() case AltHold_MotorStopped: attitude_control->reset_rate_controller_I_terms(); - attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index bc70018062..fedf1b8231 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -50,14 +50,14 @@ void ModeStabilize_Heli::run() switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: // Motors Stopped - attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_yaw_target_and_rate(false); attitude_control->reset_rate_controller_I_terms(); break; case AP_Motors::SpoolState::GROUND_IDLE: // If aircraft is landed, set target heading to current and reset the integrator // Otherwise motors could be at ground idle for practice autorotation if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) { - attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_yaw_target_and_rate(false); attitude_control->reset_rate_controller_I_terms_smoothly(); } break;