mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
eased up on the i term blocker
This commit is contained in:
parent
f71949de2e
commit
64cb2a54cf
@ -121,7 +121,8 @@ get_nav_throttle(int32_t z_error)
|
||||
{
|
||||
int16_t rate_error;
|
||||
|
||||
float dt = (abs(z_error) < 200) ? .1 : 0.0;
|
||||
float dt = (abs(z_error) < 400) ? .1 : 0.0;
|
||||
//float dt = .1;
|
||||
|
||||
// limit error to prevent I term run up
|
||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
||||
|
Loading…
Reference in New Issue
Block a user