mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
b6bd5b77c5
|
@ -187,7 +187,7 @@ get_nav_throttle(int32_t z_error)
|
|||
output = constrain((int)g.pi_throttle.get_p(rate_error), -160, 180);
|
||||
|
||||
// a positive climb rate means we're going up
|
||||
rate_d = ((rate_d + climb_rate)>>1) * 1; // replace with gain
|
||||
rate_d = ((rate_d + climb_rate)>>1) * .1; // replace with gain
|
||||
|
||||
// slight adjustment to alt hold output
|
||||
output -= constrain(rate_d, -25, 25);
|
||||
|
|
Loading…
Reference in New Issue