Upped some gains on alt hold based on testing.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3280 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-09-05 18:52:26 +00:00
parent 90187e2859
commit dd392f8c0a
1 changed files with 1 additions and 1 deletions

View File

@ -1201,7 +1201,7 @@ void update_throttle_mode(void)
case THROTTLE_AUTO:
if(invalid_throttle){
// get the AP throttle
nav_throttle = get_nav_throttle(altitude_error, 150); //150 = target speed of 1.5m/s
nav_throttle = get_nav_throttle(altitude_error, 200); //150 = target speed of 1.5m/s
// apply throttle control
g.rc_3.servo_out = get_throttle(nav_throttle);