mirror of https://github.com/ArduPilot/ardupilot
ACM: system.pde - removed reset_nav_I() to consolidate the wind control reset.
This commit is contained in:
parent
92ff8a75d5
commit
e42c64f94e
|
@ -532,8 +532,6 @@ static void set_mode(byte mode)
|
||||||
reset_nav_params();
|
reset_nav_params();
|
||||||
// remove the wind compenstaion
|
// remove the wind compenstaion
|
||||||
reset_wind_I();
|
reset_wind_I();
|
||||||
// Clears the WP navigation speed compensation
|
|
||||||
reset_nav_I();
|
|
||||||
// Clears the alt hold compensation
|
// Clears the alt hold compensation
|
||||||
reset_throttle_I();
|
reset_throttle_I();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue