diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index ba75827fca..c228f45035 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -273,18 +273,6 @@ static void throttle_slew_limit() } -// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc. -// Keeps outdated data out of our calculations -static void reset_I(void) -{ - g.pidNavRoll.reset_I(); - g.pidNavPitchAirspeed.reset_I(); - g.pidNavPitchAltitude.reset_I(); - g.pidTeThrottle.reset_I(); - g.pidWheelSteer.reset_I(); -// g.pidAltitudeThrottle.reset_I(); -} - /* We want to supress the throttle if we think we are on the ground and in an autopilot controlled throttle mode. Disable throttle if following conditions are met: diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index f1037049d0..2237a8458f 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -6,11 +6,6 @@ static void handle_process_nav_cmd() { - // reset navigation integrators - // ------------------------- - reset_I(); - - // set land_complete to false to stop us zeroing the throttle land_complete = false; diff --git a/ArduPlane/control_modes.pde b/ArduPlane/control_modes.pde index d21bc8dfdc..a8eabfa076 100644 --- a/ArduPlane/control_modes.pde +++ b/ArduPlane/control_modes.pde @@ -33,10 +33,6 @@ static void read_control_switch() oldSwitchPosition = switchPosition; prev_WP = current_loc; - - // reset navigation integrators - // ------------------------- - reset_I(); } if (g.reset_mission_chan != 0 && diff --git a/ArduPlane/events.pde b/ArduPlane/events.pde index f248fc2bd9..f863719e7c 100644 --- a/ArduPlane/events.pde +++ b/ArduPlane/events.pde @@ -75,10 +75,6 @@ static void failsafe_short_off_event() (g.short_fs_action == 1 && control_mode == RTL)) { reset_control_switch(); } - - // Reset control integrators - // --------------------- - reset_I(); } #if BATTERY_EVENT == ENABLED diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 98dcbfd6c8..cb027140f6 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -25,6 +25,12 @@ PID::get_pid(int32_t error, float scaler) if (_last_t == 0 || dt > 1000) { dt = 0; + + // if this PID hasn't been used for a full second then zero + // the intergator term. This prevents I buildup from a + // previous fight mode from causing a massive return before + // the integrator gets a chance to correct itself + _integrator = 0; } _last_t = tnow;