mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-13 03:18:29 -04:00
temp removed alt D term until more testing
This commit is contained in:
parent
e6ec80bb21
commit
f25d741f62
@ -187,10 +187,10 @@ get_nav_throttle(int32_t z_error)
|
|||||||
output = constrain((int)g.pi_throttle.get_p(rate_error), -160, 180);
|
output = constrain((int)g.pi_throttle.get_p(rate_error), -160, 180);
|
||||||
|
|
||||||
// a positive climb rate means we're going up
|
// 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
|
// slight adjustment to alt hold output
|
||||||
output -= constrain(rate_d, -25, 25);
|
//output -= constrain(rate_d, -25, 25);
|
||||||
|
|
||||||
// light filter of output
|
// light filter of output
|
||||||
output = (old_output * 3 + output) / 4;
|
output = (old_output * 3 + output) / 4;
|
||||||
|
Loading…
Reference in New Issue
Block a user