mirror of https://github.com/ArduPilot/ardupilot
made resetting throttle cruise a function
This commit is contained in:
parent
589f8bc557
commit
c970ba4f93
|
@ -1877,17 +1877,11 @@ 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.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
|
||||
update_throttle_cruise();
|
||||
}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.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
|
||||
update_throttle_cruise();
|
||||
}else {
|
||||
manual_boost = 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue