mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM: Attitude.pde - consolidated wind I term resets
This commit is contained in:
parent
e42c64f94e
commit
722a4d01e8
@ -255,7 +255,6 @@ static void reset_I_all(void)
|
||||
{
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
reset_nav_I();
|
||||
reset_wind_I();
|
||||
reset_throttle_I();
|
||||
reset_optflow_I();
|
||||
@ -282,13 +281,14 @@ static void reset_optflow_I(void)
|
||||
static void reset_wind_I(void)
|
||||
{
|
||||
// Wind Compensation
|
||||
// this i is not currently being used, but we reset it anyway
|
||||
// because someone may modify it and not realize it, causing a bug
|
||||
g.pi_loiter_lat.reset_I();
|
||||
g.pi_loiter_lon.reset_I();
|
||||
}
|
||||
|
||||
static void reset_nav_I(void)
|
||||
{
|
||||
// Rate control for WP navigation
|
||||
g.pid_loiter_rate_lat.reset_I();
|
||||
g.pid_loiter_rate_lon.reset_I();
|
||||
|
||||
g.pid_nav_lat.reset_I();
|
||||
g.pid_nav_lon.reset_I();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user