From 63f8491ad3c58f8b45e6c60453a36eb30acc0da9 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Mon, 28 Mar 2011 16:11:08 +0000 Subject: [PATCH] RC_3 - the throttle channel dead zone upped to 60 to avoid noise issues git-svn-id: https://arducopter.googlecode.com/svn/trunk@1825 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/radio.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopterMega/radio.pde b/ArduCopterMega/radio.pde index 371a69f7a1..4b837f86d1 100644 --- a/ArduCopterMega/radio.pde +++ b/ArduCopterMega/radio.pde @@ -19,7 +19,7 @@ void init_rc_in() // set rc dead zones g.rc_1.dead_zone = 60; // 60 = .6 degrees g.rc_2.dead_zone = 60; - g.rc_3.dead_zone = 20; + g.rc_3.dead_zone = 60; g.rc_4.dead_zone = 500; //set auxiliary ranges