From dd392f8c0a74fa0ff603ae5283792cd335fcdfcb Mon Sep 17 00:00:00 2001 From: jasonshort Date: Mon, 5 Sep 2011 18:52:26 +0000 Subject: [PATCH] Upped some gains on alt hold based on testing. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3280 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/ArduCopterMega.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopterMega/ArduCopterMega.pde b/ArduCopterMega/ArduCopterMega.pde index 6a4afefeb1..f89b9ffb8f 100644 --- a/ArduCopterMega/ArduCopterMega.pde +++ b/ArduCopterMega/ArduCopterMega.pde @@ -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);