mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
Alt hold fix
This commit is contained in:
parent
c7ac328613
commit
0446cae242
@ -94,12 +94,10 @@ get_nav_throttle(long z_error)
|
|||||||
// limit error to prevent I term run up
|
// limit error to prevent I term run up
|
||||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
||||||
int rate_error = g.pi_alt_hold.get_pi(z_error, .1); //_p = .85
|
int rate_error = g.pi_alt_hold.get_pi(z_error, .1); //_p = .85
|
||||||
|
|
||||||
rate_error = rate_error - climb_rate;
|
rate_error = rate_error - climb_rate;
|
||||||
|
|
||||||
// limit the rate
|
// limit the rate
|
||||||
rate_error = constrain(rate_error, -80, 140);
|
return constrain((int)g.pi_throttle.get_pi(rate_error, .1), -120, 180);
|
||||||
return (int)g.pi_throttle.get_pi(rate_error, .1);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static int
|
static int
|
||||||
|
Loading…
Reference in New Issue
Block a user