mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Altitude hold bug fix - changed g.throttle_cruise to be updated to steal I term from correct controller
This commit is contained in:
parent
156b496bab
commit
755cb4b201
@ -1280,14 +1280,14 @@ adjust_altitude()
|
||||
// we remove 0 to 100 PWM from hover
|
||||
manual_boost = g.rc_3.control_in - 180;
|
||||
manual_boost = max(-120, manual_boost);
|
||||
g.throttle_cruise += g.pi_alt_hold.get_integrator();
|
||||
g.throttle_cruise += g.pi_throttle.get_integrator();
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
|
||||
}else if (g.rc_3.control_in >= 650){
|
||||
// we add 0 to 100 PWM to hover
|
||||
manual_boost = g.rc_3.control_in - 650;
|
||||
g.throttle_cruise += g.pi_alt_hold.get_integrator();
|
||||
g.throttle_cruise += g.pi_throttle.get_integrator();
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user