From 470a60f8284aff59a462eff57179846ecf3c8f99 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 22 Aug 2019 20:07:43 +1000 Subject: [PATCH] Plane: reset steering in MANUAL or when not stabilising --- ArduPlane/Attitude.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index febda075be..465eb61da6 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -363,7 +363,9 @@ void Plane::stabilize_acro(float speed_scaler) void Plane::stabilize() { if (control_mode == &mode_manual) { - // nothing to do + // reset steering controls + steer_state.locked_course = false; + steer_state.locked_course_err = 0; return; } float speed_scaler = get_speed_scaler(); @@ -384,6 +386,10 @@ void Plane::stabilize() rollController.reset_I(); pitchController.reset_I(); yawController.reset_I(); + + // and reset steering controls + steer_state.locked_course = false; + steer_state.locked_course_err = 0; } last_stabilize_ms = now;