AltHold - another correction to the manual boost. Hopefully properly transferring building up I terms to g.throttle_cruise

This commit is contained in:
unknown 2011-11-06 19:06:13 +08:00
parent 28032d0561
commit 8ca8ca3e73

View File

@ -1284,14 +1284,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_throttle.get_integrator();
g.throttle_cruise += (g.pi_alt_hold.get_integrator() * g.pi_throttle.kP() + 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_throttle.get_integrator();
g.throttle_cruise += (g.pi_alt_hold.get_integrator() * g.pi_throttle.kP() + g.pi_throttle.get_integrator());
g.pi_alt_hold.reset_I();
g.pi_throttle.reset_I();