diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index f475e7ffc8..885772e66f 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -541,6 +541,8 @@ void Mode::make_safe_ground_handling(bool force_throttle_unlimited) break; } + pos_control->relax_velocity_controller_xy(); + pos_control->update_xy_controller(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero pos_control->update_z_controller(); // we may need to move this out diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index f3b084491f..25d6942f80 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -892,7 +892,6 @@ void ModeAuto::wp_run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - wp_nav->wp_and_spline_init(); return; } @@ -989,7 +988,6 @@ void ModeAuto::loiter_run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - wp_nav->wp_and_spline_init(); return; } @@ -1015,7 +1013,7 @@ void ModeAuto::loiter_to_alt_run() { // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately if (is_disarmed_or_landed() || !motors->get_interlock()) { - zero_throttle_and_relax_ac(); + make_safe_ground_handling(); return; } diff --git a/ArduCopter/mode_brake.cpp b/ArduCopter/mode_brake.cpp index dae8ecdb65..55d71f1c63 100644 --- a/ArduCopter/mode_brake.cpp +++ b/ArduCopter/mode_brake.cpp @@ -37,7 +37,6 @@ void ModeBrake::run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - pos_control->relax_velocity_controller_xy(); pos_control->relax_z_controller(0.0f); return; }