APM: reset steering PID integrator in reset_I()
This commit is contained in:
parent
3d0ef1b3e6
commit
9fbdcdcf84
@ -273,6 +273,7 @@ static void reset_I(void)
|
|||||||
g.pidNavPitchAirspeed.reset_I();
|
g.pidNavPitchAirspeed.reset_I();
|
||||||
g.pidNavPitchAltitude.reset_I();
|
g.pidNavPitchAltitude.reset_I();
|
||||||
g.pidTeThrottle.reset_I();
|
g.pidTeThrottle.reset_I();
|
||||||
|
g.pidWheelSteer.reset_I();
|
||||||
// g.pidAltitudeThrottle.reset_I();
|
// g.pidAltitudeThrottle.reset_I();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user