mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
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:
parent
d93861f4d2
commit
d13d117e61
@ -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.
|
/* 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:
|
Disable throttle if following conditions are met:
|
||||||
|
@ -6,11 +6,6 @@
|
|||||||
static void
|
static void
|
||||||
handle_process_nav_cmd()
|
handle_process_nav_cmd()
|
||||||
{
|
{
|
||||||
// reset navigation integrators
|
|
||||||
// -------------------------
|
|
||||||
reset_I();
|
|
||||||
|
|
||||||
|
|
||||||
// set land_complete to false to stop us zeroing the throttle
|
// set land_complete to false to stop us zeroing the throttle
|
||||||
land_complete = false;
|
land_complete = false;
|
||||||
|
|
||||||
|
@ -33,10 +33,6 @@ static void read_control_switch()
|
|||||||
|
|
||||||
oldSwitchPosition = switchPosition;
|
oldSwitchPosition = switchPosition;
|
||||||
prev_WP = current_loc;
|
prev_WP = current_loc;
|
||||||
|
|
||||||
// reset navigation integrators
|
|
||||||
// -------------------------
|
|
||||||
reset_I();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (g.reset_mission_chan != 0 &&
|
if (g.reset_mission_chan != 0 &&
|
||||||
|
@ -75,10 +75,6 @@ static void failsafe_short_off_event()
|
|||||||
(g.short_fs_action == 1 && control_mode == RTL)) {
|
(g.short_fs_action == 1 && control_mode == RTL)) {
|
||||||
reset_control_switch();
|
reset_control_switch();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Reset control integrators
|
|
||||||
// ---------------------
|
|
||||||
reset_I();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if BATTERY_EVENT == ENABLED
|
#if BATTERY_EVENT == ENABLED
|
||||||
|
@ -25,6 +25,12 @@ PID::get_pid(int32_t error, float scaler)
|
|||||||
|
|
||||||
if (_last_t == 0 || dt > 1000) {
|
if (_last_t == 0 || dt > 1000) {
|
||||||
dt = 0;
|
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;
|
_last_t = tnow;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user