More power to descend

This commit is contained in:
Jason Short 2011-12-15 16:09:44 -08:00
parent bfab9f52e9
commit 4e280bb0dc
1 changed files with 2 additions and 2 deletions

View File

@ -121,7 +121,7 @@ get_stabilize_yaw(int32_t target_angle)
return (int)rate + iterm;
}
#define ALT_ERROR_MAX 300
#define ALT_ERROR_MAX 400
static int16_t
get_nav_throttle(int32_t z_error)
{
@ -143,7 +143,7 @@ get_nav_throttle(int32_t z_error)
rate_error = rate_error - climb_rate;
// limit the rate
rate_error = constrain((int)g.pi_throttle.get_pi(rate_error, .1), -120, 180);
rate_error = constrain((int)g.pi_throttle.get_pi(rate_error, .1), -160, 180);
// output control:
return rate_error + iterm;