APM: removed reset_I() and instead auto-reset integrator in PID library

this prevents us resetting key integrators on waypoint change, while
still preventing old integrators being used when a PID starts to be
used again
This commit is contained in:
Andrew Tridgell 2012-08-27 16:58:40 +10:00
parent 93cde71180
commit fc942b2ff9
5 changed files with 6 additions and 25 deletions

View File

@ -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:

View File

@ -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;

View File

@ -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 &&

View File

@ -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

View File

@ -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;