mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
removed debugging code
This commit is contained in:
parent
d5fb801678
commit
ccc2746a22
@ -94,7 +94,7 @@ get_nav_throttle(int32_t z_error)
|
||||
bool calc_i = (abs(z_error) < ALT_ERROR_MAX);
|
||||
// limit error to prevent I term run up
|
||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
||||
int rate_error = g.pi_alt_hold.get_pi(z_error, .1, false); //_p = .85
|
||||
int rate_error = g.pi_alt_hold.get_pi(z_error, .1, calc_i); //_p = .85
|
||||
rate_error = rate_error - climb_rate;
|
||||
|
||||
// limit the rate
|
||||
|
Loading…
Reference in New Issue
Block a user