mirror of https://github.com/ArduPilot/ardupilot
ACM: increased the available rate error constrain, it was too low
This commit is contained in:
parent
285f2dd791
commit
bb56cea1ac
|
@ -192,7 +192,7 @@ get_nav_throttle(int32_t z_error)
|
|||
|
||||
// convert to desired Rate:
|
||||
rate_error = g.pi_alt_hold.get_p(z_error);
|
||||
rate_error = constrain(rate_error, -150, 150);
|
||||
rate_error = constrain(rate_error, -250, 250);
|
||||
|
||||
// limit error to prevent I term wind up
|
||||
z_error = constrain(z_error, -400, 400);
|
||||
|
|
Loading…
Reference in New Issue