mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
increased the rate error for more responsive alt hold
This commit is contained in:
parent
a924c3685e
commit
1ce267f904
@ -203,7 +203,7 @@ get_nav_throttle(int32_t z_error)
|
|||||||
|
|
||||||
// convert to desired Rate:
|
// convert to desired Rate:
|
||||||
rate_error = g.pi_alt_hold.get_p(z_error);
|
rate_error = g.pi_alt_hold.get_p(z_error);
|
||||||
rate_error = constrain(rate_error, -100, 100);
|
rate_error = constrain(rate_error, -150, 150);
|
||||||
|
|
||||||
// limit error to prevent I term wind up
|
// limit error to prevent I term wind up
|
||||||
z_error = constrain(z_error, -400, 400);
|
z_error = constrain(z_error, -400, 400);
|
||||||
|
Loading…
Reference in New Issue
Block a user