diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index 0fd6148c5a..b8c33bd657 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -56,9 +56,6 @@ bool Mode::enter() plane.auto_state.vtol_mode = false; plane.auto_state.vtol_loiter = false; - // reset steering integrator on mode change - plane.steerController.reset_I(); - bool enter_result = _enter(); if (enter_result) { @@ -69,6 +66,12 @@ bool Mode::enter() plane.throttle_suppressed = plane.auto_throttle_mode; plane.adsb.set_is_auto_mode(plane.auto_navigation_mode); + + // reset steering integrator on mode change + plane.steerController.reset_I(); + + // update RC failsafe, as mode change may have necessitated changing the failsafe throttle + plane.control_failsafe(); } return enter_result; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 304ba7ff68..b74587176f 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -260,25 +260,11 @@ bool Plane::set_mode(Mode &new_mode, const mode_reason_t reason) previous_mode_reason = control_mode_reason; control_mode_reason = reason; -#if CAMERA == ENABLED - camera.set_is_auto_mode(control_mode == &mode_auto); -#endif - if (previous_mode == &mode_autotune && control_mode != &mode_autotune) { // restore last gains autotune_restore(); } - // zero initial pitch and highest airspeed on mode change - auto_state.highest_airspeed = 0; - auto_state.initial_pitch_cd = ahrs.pitch_sensor; - - // disable taildrag takeoff on mode change - auto_state.fbwa_tdrag_takeoff_mode = false; - - // start with previous WP at current location - prev_WP_loc = current_loc; - // attempt to enter new mode if (!new_mode.enter()) { // Log error that we failed to enter desired flight mode @@ -301,12 +287,6 @@ bool Plane::set_mode(Mode &new_mode, const mode_reason_t reason) logger.Write_Mode(control_mode->mode_number(), control_mode_reason); notify_mode(*control_mode); - // reset steering integrator on mode change - steerController.reset_I(); - - // update RC failsafe, as mode change may have necessitated changing the failsafe throttle - control_failsafe(); - return true; }